Skip to content

ArduPlane: enable soaring in LOITER and GUIDED modes#32034

Open
Maarrk wants to merge 2 commits into
ArduPilot:masterfrom
Maarrk:pr-soaring-modes
Open

ArduPlane: enable soaring in LOITER and GUIDED modes#32034
Maarrk wants to merge 2 commits into
ArduPilot:masterfrom
Maarrk:pr-soaring-modes

Conversation

@Maarrk
Copy link
Copy Markdown
Contributor

@Maarrk Maarrk commented Jan 27, 2026

  • Moved soaring altitude target to a function to reuse the same logic in LOITER and GUIDED modes.
  • When soaring is interrupted with a switch, FBWB, LOITER and GUIDED maintain current altitude.

These changes are motivated by practical usage of Soaring functionality in a @FlyfocusUAV airplane. We would benefit a lot from having it available when using "click on map to fly there". I understand that changes to mode behaviour should not be enabled by default, and instead controlled with some configuration. My first choice is a new FlightOption but I'd like to hear some input on that.

The behavior was tested in SITL and works as intended. The changes compile for all targets with Tools/scripts/build_all.sh, and commit was made with Tools/gittools/git-subsystems-split.

@Maarrk Maarrk marked this pull request as ready for review February 4, 2026 14:10
Comment thread ArduPlane/mode_loiter.cpp Outdated
Comment thread ArduPlane/mode_guided.cpp Outdated
Comment thread ArduPlane/navigation.cpp Outdated
Comment thread ArduPlane/soaring.cpp Outdated
@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented Feb 5, 2026

Thank you @magicrub for the quick review, I applied the suggested changes with some explanation about soaring_was_active

@Maarrk Maarrk requested a review from magicrub February 5, 2026 11:24
@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Feb 5, 2026
@IamPete1
Copy link
Copy Markdown
Member

Its not clear why the goal is here, you explain very well what the PR does but not the why, what is the extra functionality that this change gives?

@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented Feb 12, 2026

We found that in practice we control the fixed-wing mostly by "click on map to fly there". Currently that is Guided mode. Endurance would improve if soaring were available there, even climb and glide without getting thermals seems to be beneficial on our glider. If there is another way to get that result, I'm happy to rework this feature, possibly with some adjustments in ground control software, but for now that's what we found.

Auto mode isn't a good solution for us, because for fixed-wing (where soaring is applicable), there is some considerable effort in planning the landing, so the operator doesn't modify the mission ad hoc.

@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented Feb 12, 2026

Re: @IamPete1 I don't think accepting target position in Thermal mode would be the same, because when there's no lift to be found the autopilot will exit this mode, and we're interested in gliding along a route as well.

Copy link
Copy Markdown
Contributor

@Georacer Georacer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The motivation of this PR and the way it's done seams reasonable to me.
I'm speaking as a non-soaring expert here, of course.

But we definitely need some new autotests for this functionality, or edits in the existing autotest for soaring.

Comment thread ArduPlane/mode_guided.cpp
#endif // AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
{
#if HAL_SOARING_ENABLED
plane.set_soaring_altitude();
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm a bit hesitant with this. In FBWB and CRUISE the pilot files VLOS or at least VLOS.
But with LOITER and GUIDED, terrain becomes an issue. How will this play nice with a terrain where ALT_CUTOFF+10+<home_alt> is still lower than the terrain elevation?

Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Perhaps an answer to my question would be "the same way this is treated in AUTO".

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

All altitudes SOAR_ALT_MIN, SOAR_ALT_CUTOFF and SOAR_ALT_MAX are relative to home. Currently there no exceptions to that, including AUTO mode.


If we were to support a terrain height check, I think we should make it follow the present Terrain Following feature. Add another bit to TERRAIN_FOLLOW for Soaring and then check SOAR_ALT_MIN against terrain instead of home if that bit is set. But I think that both regarding code and user experience that is a separate feature that we can discuss in a separate Issue/PR if you think it's a requirement for GUIDED

Copy link
Copy Markdown
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Needs an autotest

Comment thread ArduPlane/mode.h Outdated
const char *name() const override { return "Loiter"; }
const char *name4() const override { return "LOIT"; }

bool does_automatic_thermal_switch() const override { return true; }
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Move this down to the other does method declarations - similarly in other file

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There were more modes with that ordering in the same file, I moved them around as you suggested. I don't know what other file you were referring to, I'd like you to confirm this

Comment thread ArduPlane/mode_guided.cpp Outdated
Comment thread ArduPlane/mode_loiter.cpp
plane.update_fbwb_speed_height();
} else {
plane.calc_nav_pitch();
#if HAL_SOARING_ENABLED
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Copy/paste problem - make a method in the base class

Copy link
Copy Markdown
Contributor Author

@Maarrk Maarrk Feb 23, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I moved as much logic as I can to the set_soaring_altitude function of Plane, but the modes manage their internal state a bit differently, I don't think I can factor it out anymore.

Now the function has considerably more complicated return value, but it's documented at declaration and all call sites.

Comment thread ArduPlane/soaring.cpp Outdated
Comment thread ArduPlane/soaring.cpp Outdated
@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented Feb 23, 2026

@Georacer, @peterbarker I extended the existing Soaring autotest. In the section without thermals, I added the following changes related to this PR:

  • GUIDED glides and climbs when soaring is enabled
  • LOITER glides and climbs when soaring is enabled
  • All tested modes maintain current altitude when soaring is interrupted with the switch (altitude ±5m after 10s)

Verified that it succeeds on my machine with: Tools/autotest/autotest.py build.Plane test.Plane.Soaring

@Maarrk Maarrk force-pushed the pr-soaring-modes branch 2 times, most recently from 88b99bc to bed74a2 Compare February 23, 2026 09:13
@Georacer
Copy link
Copy Markdown
Contributor

@Maarrk the soaring test does seem to fail. Perhaps something slipped through?

…de on exit.

Co-authored-by: Julian <53869112+zyromskij@users.noreply.github.com>
Reviewed-by: Peter Barker <pbarker@barker.dropbear.id.au>
@Maarrk Maarrk force-pushed the pr-soaring-modes branch from bed74a2 to 6bb4edd Compare March 2, 2026 09:38
…n exit.

Co-authored-by: Julian <53869112+zyromskij@users.noreply.github.com>
Reviewed-by: Peter Barker <pbarker@barker.dropbear.id.au>
@Maarrk Maarrk force-pushed the pr-soaring-modes branch from 6bb4edd to a77258e Compare March 2, 2026 09:46
@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented Mar 2, 2026

It turns out that the simulation hit terrain at 62m relative altitude. Probably an unfortunate timing of exiting some circling towards a mountain. I fixed it by increasing SOAR_ALT_MIN above that height (which a regular user should do in mountainous terrain).

Also adjusted the "maintain altitude when disabling soaring" checks to wait longer but have a wider altitude tolerance, for more repeatable tests.

Copy link
Copy Markdown
Contributor

@Georacer Georacer left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this PR indeed does what it advertises and doesn't break existing functionality.

BUT it really needs the corresponding wiki changes. The introduced functionality, albeit useful is a bit complex and needs good documentation.

Comment thread ArduPlane/navigation.cpp
// Just stopped soaring in this mode

// Continue flying with current altitude
plane.set_target_altitude_current();
Copy link
Copy Markdown
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let me see if I get this right.

Before:

  • If soaring was active
    • and throttle was suppressed, we would maintain altitude.
    • otherwise we would climb to min soaring alt.
  • Otherwise do nothing.

Now:

  • (entering set_soaring_altitude()) If soaring is not active, then return True the first time.
    • Set the altitude target to the current altitude.
    • The second time over, nothing will happen. Alt. control goes as usual.
  • If soaring is active
    • and throttle is suppressed, then let altitude glide down.
    • otherwise climb to min soaring alt.
    • FINALLY return false (returned to update_fbwb_speed_height() and do nothing more.

It's a bit complicated, but right now I don't have an alternative at hand.

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Before:

If soaring was active
and throttle was suppressed, we would maintain altitude.

We would actually let the aircraft glide down, since throttle is suppressed.

otherwise we would climb to min soaring alt.

This code was moved to set_soaring_altitude because previously the same logic was in a bunch of places.

I know this call site got a bit more involved, but on the request of @peterbarker now the switching logic is provided from only one place. The return value of the function is there to allow the mode calling it to know "we just ended soaring". I couldn't do the "maintain current altitude" feature from soaring itself, because it's a bit different for each supported flight mode. Most importantly, the behaviour is not complicated from end user's perspective:

In supported modes (not AUTO) the vehicle will maintain current altitude when soaring is disabled.
quoted from ArduPilot/ardupilot_wiki#7457)

I feel that this is easy to understand, but also makes sense that we don't lose all the energy we saved on powered climb to what FBWB happened to be flying before a thermal was detected.


BUT it really needs the corresponding wiki changes.

Completely agree, and I think it would be fair to introduce "Merge on wiki completion" policy for user-facing features. But that's a discussion for another day :)

@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented May 6, 2026

The wiki is written in ArduPilot/ardupilot_wiki#7457, I believe I already addressed all code suggestions, can I get some update what's blocking the merge?

@rmackay9
Copy link
Copy Markdown
Contributor

rmackay9 commented May 6, 2026

Hi @Maarrk, I've added it to the DevCall agenda so it'll at least be reviewed then

@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented May 8, 2026

@rmackay9 if you mean the call on 2026-05-11, that starts on my midnight but I'll see if I manage to attend. Thanks for your consideration!

@rmackay9
Copy link
Copy Markdown
Contributor

rmackay9 commented May 8, 2026

Hi @Maarrk,

Alternatively we could add it to the EUDevCall which is at 4pm JST time on Wednesdays. The timing of the dev calls is on this wiki page.

@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented May 9, 2026

Thanks @rmackay9, but funnily enough Wednesday morning doesn't work for me, I'll see you on Monday with caffeine by my side

Copy link
Copy Markdown
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we should add a soaring parameter with bits (maybe even the enable param) to enable/disable soaring in these modes. If I understand correctly once this is merged everyone with soaring enabled will get soaring in loiter and guided if they want it or not.

Comment thread ArduPlane/mode_loiter.cpp
Comment on lines +37 to +38
plane.set_target_altitude_current();
plane.next_WP_loc.set_alt_cm(plane.target_altitude.amsl_cm, Location::AltFrame::ABSOLUTE);
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't think this will work correctly if terrain following is enabled? I see we follow the same pattern for nav-scripting, but that might well be wrong too.

To test make sure that terrain following works before and after soaring kicks in.

Copy link
Copy Markdown
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I haven't done any work with terrain following, I will familiarise myself with this feature and test/autotest it, thanks for the hint

Comment thread ArduPlane/soaring.cpp
// through SOAR_ALT_CUTOFF, thus triggering throttle suppression and return to glide.
target_altitude.amsl_cm = 100 * (plane.g2.soaring_controller.get_alt_cutoff() + 10) + AP::ahrs().get_home().alt;
}
soaring_was_active = true;
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This flag is only kept upto date in the new modes, it needs to be cleared when changing to a mode that does not support soaring. Maybe clear it in the init_cruising function?

@Maarrk
Copy link
Copy Markdown
Contributor Author

Maarrk commented May 11, 2026

I think we should add a soaring parameter with bits (maybe even the enable param) to enable/disable soaring in these modes. If I understand correctly once this is merged everyone with soaring enabled will get soaring in loiter and guided if they want it or not.

Your understanding is correct @IamPete1, I agree we should put it behind some bitmask:

I understand that changes to mode behaviour should not be enabled by default, and instead controlled with some configuration. My first choice is a new FlightOption but I'd like to hear some input on that.

@rmackay9
Copy link
Copy Markdown
Contributor

Hi @Maarrk, we briefly discussed this at the dev call but we decided you already had some feedback from @IamPete1 to take care of. Feel free to ping us again if it gets stuck and we can add it back to the call

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

WikiNeeded needs wiki update

Projects

Status: No status

Development

Successfully merging this pull request may close these issues.

8 participants